39d9520edd48a02f8dac2ebda117529bddad065c,TeamCode/src/main/java/org/firstinspires/ftc/teamcode/JellyfishTeleopOmni_Linear.java,JellyfishTeleopOmni_Linear,runOpMode,#,45
Before Change
}
if (gamepad2.dpad_up && gamepad2.left_trigger > 0) {
leftflywheelSpeed -= FLYWHEEL_SPEED_INCREMENT;
leftflywheelSpeed = Range.clip(leftflywheelSpeed, INITIAL_FLYWHEEL_SPEED, 1.0);
robot.flywheelLeftMotorRampControl.setPowerTo(leftflywheelSpeed);
//
// }
//motors start slow and get faster
robot.flywheelLeftMotorRampControl.checkMotor();
robot.flywheelRightMotorRampControl.checkMotor();
// Send telemetry message to signify robot running;
telemetry.addData("Clear", robot.colorSensor.alpha());
telemetry.addData("Red ", robot.colorSensor.red());
telemetry.addData("Green", robot.colorSensor.green());
telemetry.addData("Blue ", robot.colorSensor.blue());
telemetry.addData("Raw Left", "%.2f", robot.odsSensorL.getRawLightDetected());
telemetry.addData("Raw Right", "%.2f", robot.odsSensorR.getRawLightDetected());
telemetry.addData("Y", "%.2f", gamepad1.right_stick_y);
telemetry.addData("X", "%.2f", gamepad1.right_stick_x);
//telemetry.addData("Hue", hsvValues[0]);
//telemetry.addData("conveyer", "%.2f", robot.conveyerBeltMotor.getPower());
telemetry.addData("gyro", "%7d", robot.gyro.getHeading());
telemetry.update();
After Change
}
if (gamepad2.dpad_up && gamepad2.left_bumper) {
leftflywheelSpeed -= FLYWHEEL_SPEED_INCREMENT;
leftflywheelSpeed = Range.clip(leftflywheelSpeed, INITIAL_FLYWHEEL_SPEED, 1.0);
robot.flywheelLeftMotorRampControl.setPowerTo(leftflywheelSpeed);
}
//motors start slow and get faster
robot.flywheelLeftMotorRampControl.checkMotor();
// robot.flywheelRightMotorRampControl.checkMotor();
// Send telemetry message to signify robot running;
telemetry.addData("Clear", robot.colorSensor.alpha());
telemetry.addData("Red ", robot.colorSensor.red());
telemetry.addData("Green", robot.colorSensor.green());
telemetry.addData("Blue ", robot.colorSensor.blue());
telemetry.addData("Raw Left", "%.2f", robot.odsSensorL.getRawLightDetected());
telemetry.addData("Raw Right", "%.2f", robot.odsSensorR.getRawLightDetected());
telemetry.addData("Y", "%.2f", gamepad1.right_stick_y);
telemetry.addData("X", "%.2f", gamepad1.right_stick_x);
//telemetry.addData("Hue", hsvValues[0]);
telemetry.addData("gyro", "%7d", robot.gyro.getHeading());
telemetry.update();